7. Rigorous error bounds using IntervalArithmetic

This example is also available as a Jupyter notebook that can be run locally The notebook can be found in the examples directory of the package. If the notebooks are missing, you may need to run using Pkg; Pkg.build().

Floating-point error

In computers, real numbers are commonly approximated using floating-point numbers, such as Julia's Float64. Unfortunately, not all real numbers can be exactly represented as a finite-size floating-point number, and the results of operations on floating-point numbers can only approximate the results of applying the operation to a true real number. This results in peculiarities like:

2.6 - 0.7 - 1.9
2.220446049250313e-16

IntervalArithmetic.jl can be used to quantify floating point error, by computing rigorous worst-case bounds on floating point error, within which the true result is guaranteed to lie.

using IntervalArithmetic
 Activating environment at `~/work/RigidBodyDynamics.jl/RigidBodyDynamics.jl/examples/7. Rigorous error bounds using IntervalArithmetic/Project.toml`

IntervalArithmetic.jl provides the Interval type, which stores an upper and a lower bound:

i = Interval(1.0, 2.0)
[1, 2]
dump(i)
IntervalArithmetic.Interval{Float64}
  lo: Float64 1.0
  hi: Float64 2.0

IntervalArithmetic.jl provides overloads for most common Julia functions that take these bounds into account. For example:

i + i
[2, 4]
sin(i)
[0.84147, 1]

Note that the bounds computed by IntervalArithmetic.jl take floating point error into account. Also note that a given real number, once converted to (approximated by) a floating-point number may not be equal to the original real number. To rigorously construct an Interval that contains a given real number as an input, IntervalArithmetic.jl provides the @interval macro:

i = @interval(2.9)
i.lo === i.hi
false
dump(i)
IntervalArithmetic.Interval{Float64}
  lo: Float64 2.9
  hi: Float64 2.9000000000000004

Compare this to

i = Interval(2.9)
i.lo === i.hi
true
dump(i)
IntervalArithmetic.Interval{Float64}
  lo: Float64 2.9
  hi: Float64 2.9

As an example, consider again the peculiar result from before, now using interval arithmetic:

i = @interval(2.6) - @interval(0.7) - @interval(1.9)
[-6.66134e-16, 2.22045e-16]

showing that the true result, 0, is indeed in the guaranteed interval, and indeed:

using Test
@test (2.6 - 0.7 - 1.9) ∈ i
Test Passed

Accuracy of RigidBodyDynamics.jl's mass_matrix

Let's use IntervalArithmetic.jl to establish rigorous bounds on the accuracy of the accuracy of the mass_matrix algorithm for the Acrobot (double pendulum) in a certain configuration. Let's get started.

using RigidBodyDynamics

We'll create a Mechanism by parsing the Acrobot URDF, passing in Interval{Float64} as the type used to store the parameters (inertias, link lengths, etc.) of the mechanism. Note that the parameters parsed from the URDF are treated as floating point numbers (i.e., like Interval(2.9) instead of @interval(2.9) above).

const T = Interval{Float64}
srcdir = dirname(pathof(RigidBodyDynamics))
urdf = joinpath(srcdir, "..", "test", "urdf", "Acrobot.urdf")
const mechanism = parse_urdf(urdf; scalar_type=T)
state = MechanismState(mechanism)
MechanismState{IntervalArithmetic.Interval{Float64}, IntervalArithmetic.Interval{Float64}, IntervalArithmetic.Interval{Float64}, …}(…)

Let's set the initial joint angle of the shoulder joint to the smallest Interval{Float64} containing the real number $1$, and similarly for the elbow joint:

shoulder, elbow = joints(mechanism)
set_configuration!(state, shoulder, @interval(1))
set_configuration!(state, elbow, @interval(2));

And now we can compute the mass matrix as normal:

M = mass_matrix(state)
2×2 LinearAlgebra.Symmetric{IntervalArithmetic.Interval{Float64},Array{IntervalArithmetic.Interval{Float64},2}}:
 [1.8307, 1.83071]     [0.913853, 0.913854]
 [0.913853, 0.913854]  [1.32999, 1.33001]

Woah, those bounds look pretty big. RigidBodyDynamics.jl must not be very accurate! Actually, things aren't so bad; the issue is just that IntervalArithmetic.jl isn't kidding when it comes to guaranteed bounds, and that includes printing the numbers in shortened form. Here are the lengths of the intervals:

err = map(x -> x.hi - x.lo, M)
2×2 Array{Float64,2}:
 3.9968e-15   4.88498e-15
 4.88498e-15  6.43929e-15
@test maximum(abs, err) ≈ 0 atol = 1e-14
Test Passed

Rigorous (worst-case) uncertainty propagation

IntervalArithmetic.jl can also be applied to propagate uncertainty in a rigorous way when the inputs themselves are uncertain. Consider for example the case that we only know the joint angles up to $\pm 0.05$ radians:

set_configuration!(state, shoulder, @interval(0.95, 1.05))
set_configuration!(state, elbow, @interval(1.95, 2.05));

and let's compute bounds on the center of mass position:

center_of_mass(state)
Point3D in "world": IntervalArithmetic.Interval{Float64}[[-0.770193, -0.630851], [0.199999, 0.200001], [0.0167304, 0.163822]]

Note that the bounds on the $y$-coordinate are very tight, since our mechanism only lives in the $x$-$z$ plane.


This page was generated using Literate.jl.